Change MAVLink function mask back to 256 (#489)
[betaflight.git] / docs / Board - CC3D.md
blobd96abce5e1f17069a5547b2465fd474534b38cb4
1 # Board - CC3D
3 The OpenPilot Copter Control 3D aka CC3D is a board more tuned to Acrobatic flying or GPS based
4 auto-piloting.  It only has one sensor, the MPU6000 SPI based Accelerometer/Gyro.
5 It also features a 16Mbit SPI based EEPROM chip.  It has 6 ports labeled as inputs (one pin each)
6 and 6 ports labeled as motor/servo outputs (3 pins each).
8 If issues are found with this board please report via the [github issue tracker](https://github.com/cleanflight/cleanflight/issues).
10 The board has a USB port directly connected to the processor.  Other boards like the Naze and Flip32
11 have an on-board USB to uart adapter which connect to the processor's serial port instead.
13 The board cannot currently be used for hexacopters/octocopters.
15 Tricopter & Airplane support is untested, please report success or failure if you try it.
17 # Pinouts
19 The 8 pin RC_Input connector has the following pinouts when used in RX_PPM/RX_SERIAL mode
21 | Pin | Function  | Notes                            |
22 | --- | --------- | -------------------------------- |
23 | 1   | Ground    |                                  |
24 | 2   | +5V       |                                  |
25 | 3   | Unused    |                                  |
26 | 4   | SoftSerial1 TX / Sonar trigger | |
27 | 5   | SoftSerial1 RX / Sonar Echo / RSSI\_ADC    | Used either for SOFTSERIAL, SONAR or RSSI\_ADC*. Only one feature can be enabled at any time. |
28 | 6   | Current   | Enable `feature CURRENT_METER`.  Connect to the output of a current sensor, 0v-3.3v input |
29 | 7   | Battery Voltage sensor | Enable `feature VBAT`. Connect to main battery using a voltage divider, 0v-3.3v input |
30 | 8   | PPM Input | Enable `feature RX_PPM` |
32 *Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input.
34 NOTE: for the CC3D\_PPM1 build PPM input is on Pin 3 and RSSI\_ADC is on Pin 8
36 The 6 pin RC_Output connector has the following pinouts when used in RX_PPM/RX_SERIAL mode
38 | Pin | Function  | Notes |
39 | --- | ----------| ------|
40 | 1   | MOTOR 1   |       |
41 | 2   | MOTOR 2   |       |
42 | 3   | MOTOR 3   |       |
43 | 4   | MOTOR 4   |       |
44 | 5   | LED Strip |       |
45 | 6   | Unused    |       |
47 The 8 pin RC_Input connector has the following pinouts when used in RX_PARALLEL_PWM mode
49 | Pin | Function | Notes |
50 | --- | ---------| ------|
51 | 1   | Ground   |       |
52 | 2   | +5V      |       |
53 | 3   | Unused   |       |
54 | 4   | CH1      |       |
55 | 5   | CH2      |       |
56 | 6   | CH3      |       |
57 | 7   | CH4/Battery Voltage sensor      | CH4 if battery voltage sensor is disabled |
58 | 8   | CH5/CH4  | CH4 if battery voltage monitor is enabled|
60 The 6 pin RC_Output connector has the following pinouts when used in RX_PARALLEL_PWM mode
62 | Pin | Function | Notes |
63 | --- | ---------| ------|
64 | 1   | MOTOR 1  |       |
65 | 2   | MOTOR 2  |       |
66 | 3   | MOTOR 3  |       |
67 | 4   | MOTOR 4  |       |
68 | 5   | Unused   |       |
69 | 6   | Unused   |       |
71 # Serial Ports
73 | Value | Identifier   | Board Markings | Notes                                     |
74 | ----- | ------------ | -------------- | ------------------------------------------|
75 | 1     | VCP          | USB PORT       |                                           |
76 | 2     | USART1       | MAIN PORT      | Connected to an MCU controllable inverter |
77 | 3     | USART3       | FLEX PORT      |                                           |
78 | 4     | SoftSerial   | RC connector   | Pins 4 and 5 (Tx and Rx respectively)     |
80 The SoftSerial port is not available when RX_PARALLEL_PWM is used. The transmission data rate is limited to 19200 baud.
82 To connect the GUI to the flight controller you just need a USB cable to use the Virtual Com Port (VCP) or you can use UART1 (Main Port).
84 CLI access is only available via the VCP by default.
86 # Main Port
88 The main port has MSP support enabled on it by default.
90 The main port is connected to an inverter which is automatically enabled as required.  For example, if the main port is used for SBus Serial RX then an external inverter is not required.
92 # Flex Port
94 The flex port will be enabled in I2C mode unless USART3 is used.  You can connect external I2C sensors and displays to this port.
96 You cannot use USART3 and I2C at the same time.
98 ## Flex port pinout
100 | Pin | Signal             | Notes                   |
101 | --- | ------------------ | ----------------------- |
102 | 1   | GND                |                         |
103 | 2   | VCC unregulated    |                         |
104 | 3   | I2C SCL / UART3 TX | 3.3v level              |
105 | 4   | I2C SDA / UART3 RX | 3.3v level (5v tolerant |
108 # Flashing
110 There are two primary ways to get INAV onto a CC3D board.
112 * Single binary image mode - best mode if you don't want to use OpenPilot.
113 * OpenPilot Bootloader compatible image mode - best mode if you want to switch between OpenPilot and INAV.
115 ## Single binary image mode.
117 The entire flash ram on the target processor is flashed with a single image.
119 The image can be flashed by using a USB to UART adapter connected to the main port when the CC3D is put into the STM32 bootloader mode, achieved by powering on the CC3D with the SBL/3.3v pads bridged.  
121 ## OpenPilot Bootloader compatible image mode.
123 The initial section of flash ram on the target process is flashed with a bootloader which can then run the code in the
124 remaining area of flash ram.
126 The OpenPilot bootloader code also allows the remaining section of flash to be reconfigured and re-flashed by the
127 OpenPilot Ground Station (GCS) via USB without requiring a USB to uart adapter.
129 The following features are not available:
130  * Display
131  * Sonar
133 # Restoring OpenPilot bootloader
135 If you have a JLink debugger, you can use JLinkExe to flash the open pilot bootloader.
137 1. Run JLinkExe `/Applications/SEGGER/JLink/JLinkExe`
138 2. `device STM32F103CB`
139 3. `r`
140 4. `h`
141 5. `loadbin opbl.bin, 0x08000000`
142 6. `q`
143 7. Re-plug CC3D.
145 Here's an example session:
148 $ /Applications/SEGGER/JLink/JLinkExe
149 SEGGER J-Link Commander V4.90c ('?' for help)
150 Compiled Aug 29 2014 09:52:38
151 DLL version V4.90c, compiled Aug 29 2014 09:52:33
152 Firmware: J-Link ARM-OB STM32 compiled Aug 22 2012 19:52:04
153 Hardware: V7.00
154 S/N: -1
155 Feature(s): RDI,FlashDL,FlashBP,JFlash,GDBFull
156 VTarget = 3.300V
157 Info: Could not measure total IR len. TDO is constant high.
158 Info: Could not measure total IR len. TDO is constant high.
159 No devices found on JTAG chain. Trying to find device on SWD.
160 Info: Found SWD-DP with ID 0x1BA01477
161 Info: Found Cortex-M3 r1p1, Little endian.
162 Info: FPUnit: 6 code (BP) slots and 2 literal slots
163 Info: TPIU fitted.
164 Cortex-M3 identified.
165 Target interface speed: 100 kHz
166 J-Link>device STM32F103CB
167 Info: Device "STM32F103CB" selected (128 KB flash, 20 KB RAM).
168 Reconnecting to target...
169 Info: Found SWD-DP with ID 0x1BA01477
170 Info: Found SWD-DP with ID 0x1BA01477
171 Info: Found Cortex-M3 r1p1, Little endian.
172 Info: FPUnit: 6 code (BP) slots and 2 literal slots
173 Info: TPIU fitted.
174 J-Link>r
175 Reset delay: 0 ms
176 Reset type NORMAL: Resets core & peripherals via SYSRESETREQ & VECTRESET bit.
177 J-Link>h
178 PC = 0800010C, CycleCnt = 00000000
179 R0 = 0000000C, R1 = 0000003F, R2 = 00000000, R3 = 00000008
180 R4 = 00003000, R5 = 023ACEFC, R6 = 200000F0, R7 = 20000304
181 R8 = 023B92BC, R9 = 00000000, R10= ED691105, R11= F626177C
182 R12= 000F0000
183 SP(R13)= 20000934, MSP= 20000934, PSP= 20000934, R14(LR) = FFFFFFFF
184 XPSR = 01000000: APSR = nzcvq, EPSR = 01000000, IPSR = 000 (NoException)
185 CFBP = 00000000, CONTROL = 00, FAULTMASK = 00, BASEPRI = 00, PRIMASK = 00
186 J-Link>loadbin opbl.bin, 0x08000000
187 Downloading file [opbl.bin]...
188 WARNING: CPU is running at low speed (8004 kHz).
189 Info: J-Link: Flash download: Flash download into internal flash skipped. Flash contents already match
190 Info: J-Link: Flash download: Total time needed: 0.898s (Prepare: 0.709s, Compare: 0.128s, Erase: 0.000s, Program: 0.000s, Verify: 0.000s, Restore: 0.059s)
191 O.K.
192 J-Link>q